Note: This tutorial assumes that you have completed the previous tutorials: Blink.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Using Time and TF

Description: This tutorial shows how to use ros::Time and TF to create a tf publisher on the Arduino.

Tutorial Level: INTERMEDIATE

Next Tutorial: Push Button

ArduinoでTFとTimeを使う

rosserial_arduinoパッケージは、roscoreのインスタンスが走っているPCやタブレットとシンクロしているArduino上でのタイムスタンプを生成するライブラリを含んでいます。このチュートリアルでは、時間にどのようにアクセスして、tfトランスフォームをパブリッシュする例を使ってみたいと思います。

コード

ArduinoのIDEのSetupのチュートリアルに従っていれば、ArduinoのIDEのメニューのros_lib->Blinkを選ぶことによって以下のスケッチを開けるはずです。

これで、以下のコードをIDEで開くはずです。

   1 /* 
   2  * rosserial Time and TF Example
   3  * Publishes a transform at current time
   4  */
   5 
   6 #include <ros.h>
   7 #include <ros/time.h>
   8 #include <tf/transform_broadcaster.h>
   9 
  10 ros::NodeHandle  nh;
  11 
  12 geometry_msgs::TransformStamped t;
  13 tf::TransformBroadcaster broadcaster;
  14 
  15 char base_link[] = "/base_link";
  16 char odom[] = "/odom";
  17 
  18 void setup()
  19 {
  20   nh.initNode();
  21   broadcaster.init(nh);
  22 }
  23 
  24 void loop()
  25 {  
  26   t.header.frame_id = odom;
  27   t.child_frame_id = base_link;
  28   t.transform.translation.x = 1.0; 
  29   t.transform.rotation.x = 0.0;
  30   t.transform.rotation.y = 0.0; 
  31   t.transform.rotation.z = 0.0; 
  32   t.transform.rotation.w = 1.0;  
  33   t.header.stamp = nh.now();
  34   broadcaster.sendTransform(t);
  35   nh.spinOnce();
  36   delay(10);
  37 }

The Code Explained

コード解説

では、コードを読み解いていきましょう。

   6 #include <ros.h>
   7 #include <ros/time.h>
   8 #include <tf/transform_broadcaster.h>
   9 

トランスフォームブロードキャスターとともに、典型的なROSの必要なものをインクルードします。

  12 geometry_msgs::TransformStamped t;
  13 tf::TransformBroadcaster broadcaster;
  14 
  15 char base_link[] = "/base_link";
  16 char odom[] = "/odom";

次に、使用するTransformStampedのメッセージとブロードキャスターをインスタンス化します。トランスフォーマーをパブリッシュする際のフレーム名を決める必要もあります。

  21   broadcaster.init(nh);

setup関数の中で、TransformBroadcasterのinit()をnodeハンドラをパラメータとして呼び出さなくてはなりません。これをしないと、ブロードキャスターが正常にパブリッシュしません。

  26   t.header.frame_id = odom;
  27   t.child_frame_id = base_link;
  28   t.transform.translation.x = 1.0; 
  29   t.transform.rotation.x = 0.0;
  30   t.transform.rotation.y = 0.0; 
  31   t.transform.rotation.z = 0.0; 
  32   t.transform.rotation.w = 1.0;  

loop関数の中で、トランスフォームのフィールド引数を埋めます。フレームIDは正しい名前にセットされて、正しい移動と回転の値がセットされます。

  33   t.header.stamp = nh.now();

nh.now()を呼ぶと、roscpp's ros::Time::now()を使ったときのように、ros::Time::now()のインスタンスとして現在の時間を返り値にします。

  34   broadcaster.sendTransform(t);
  35   nh.spinOnce();
  36   delay(10);
  37 }

最後に、トランスフォームをパブリッシュして、spinOnceを行い、またそれらを繰り返す前に少し待ちます。トランスフォームは、実際のデータからデータのフィールド変数が常に埋められますが、いつも同じ間隔でパブリッシュされるべきです。

コードを書き込む

Arduinoにコードを書き込むには、IDEの書き込み機能を使ってください。これは、他のスケッチを書き込むのと何も変わりません。

コードを実行する

さてroscoreを新しいターミナルで立ち上げてください。

roscore

次に、残りのROSにArduinoのメッセージを送り出すrosserialのクライアントアプリケーションを実行してください。正しいシリアルポートを使っているか確認してください。

rosrun rosserial_python serial_node.py /dev/ttyUSB0

最後に、トランスフォームを以下を打つことで確認できます。

rosrun tf tf_echo odom base_link

または、以下を実行しても同じです。

rosrun tf view_frames

さらに知りたいときは

Timeのインスタンスについてより詳しい情報を見るには、rosserial/Overviewをご覧ください。

Wiki: ja/rosserial_arduino/jaTutorials/Time and TF (last edited 2012-12-24 09:22:28 by Yuto Inagaki)